Note: このチュートリアルは create your own urdf file を読み終えたことを想定しています..
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using the robot state publisher on your own robot

Description: このチュートリアルでは robot state publisher を使うことで,どのようにしてロボットの状態を tf に publish できるのかを学びます.

Tutorial Level: BEGINNER

Next Tutorial: urdf と組み合わせて robot_state_publisher を使う詳しい方法は このチュートリアルを見てください

多くの関連し合う座標系を持ったロボットを扱う際に,すべてを tf に publish することは大変な作業になります.robot state publisher はこの作業を代わりにやってくれるツールです.

frames2.png

robot state publisher はロボットの状態を tf transform library に broadcast するのに役立ちます. robot state publisher は内部にロボットの運動学モデルを持っており,ロボットの Joint の位置を教えてれば robot state publisher はロボットの各 Link の3次元における位置を計算して broadcast することができます.

robot state publisher は孤立した ROS ノードとしても使えますし,ライブラリとしても使えます.

Running as a ROS node

state_publisher

robot state publisher を走らせる一番簡単な方法はノードとして使う方法です.一般ユーザにはこの方法が推奨されています. robot state publisher を走らせるには次の2つが必要です:

state_publisher のパラメータとトピックをどのように設定するかは以下のセクションをご覧ください.

Subscribed topics

joint_states (sensor_msgs/JointState)

  • joint position information

Parameters

robot_description (urdf map)

tf_prefix (string)

  • Set the tf prefix for namespace-aware publishing of transforms. See tf_prefix for more details.

publish_frequency (double)

  • Publish frequency of state publisher, default: 50Hz.

ignore_timestamp (bool)

  • If true, ignore the publish_frequency and the timestamp of joint_states and publish a tf for each of the received joint_states. Default is "false".

use_tf_static (bool)

  • Set whether to use the /tf_static latched static transform broadcaster. Default: false.

use_tf_static (bool)

  • Set whether to use the /tf_static latched static transform broadcaster. Default: true.

Example launch file

ロボットを記述した XML ファイルと Joint の位置情報のソースを設定し終えたら,次のような launch ファイルを作成してみて下さい:

  <launch>
    <node pkg="robot_state_publisher" type="state_publisher" name="rob_st_pub" >
      <remap from="robot_description" to="different_robot_description" />
      <remap from="joint_states" to="different_joint_states" />
    </node>
  </launch>

Running as a library

上級者は自作の C++ のコードからライブラリとして robot state publisher を走らせることができます.次のヘッダを include して:

  #include <robot_state_publisher/robot_state_publisher.h>

KDL tree を引数にしたコンストラクタが必要です

  RobotStatePublisher(const KDL::Tree& tree);

そして,ロボットの状態を publish したいときは毎回 publishTransforms 関数を呼んで下さい:

  // publish moving joints
  void publishTransforms(const std::map<std::string, double>& joint_positions,
                         const ros::Time& time);

  // publish fixed joints
  void publishFixedTransforms();

第一引数は Joint の名前と位置を持った map です.第二引数は Joint の位置が記録された時間です. map がすべての Joint 名を持っていなくても大丈夫です.また, 運動学モデルにはない Joint 名を持っていても構いません.しかし,運動学モデルに含まれる Joint 名を一部でも joint state publisher に伝えていないと, tf の木構造は完成しません.

Wiki: ja/robot_state_publisher/Tutorials/Using the robot state publisher on your own robot (last edited 2013-04-30 03:56:34 by EisokuKuroiwa)